A 6-axis Robotic Arm

Can engineering students turn classroom theory into real-world robotics solutions?  During my exchange program, I embarked on a journey to answer this question by building a 6-degree-of-freedom (6DOF) robotic arm.

Overview:

During my undergraduate studies in Mechanical Engineering, I undertook an exchange program in my seventh semester that offered a unique opportunity to merge academic theory with practical application. As part of this program, I designed and developed a 6DOF robotic arm -a multidisciplinary project- that integrated mechanical design, motion planning, and real-time control. Leveraging advanced tools such as ROS2 for robot communication, MoveIt2 for motion planning, and 3D printing for prototyping, I created a functional robotic system capable of precise, versatile movements. This article outlines the project’s lifecycle, from conceptualization to implementation, highlighting the engineering challenges faced and the innovative solutions employed.

Project Objectives

  1.  
    1. Gain hands-on experience with ROS2 to understand its capabilities in robot communication, control, and integration with motion planning systems.

    2. Apply forward and inverse kinematics principles to design and control the robotic arm, enhancing my knowledge of robotic motion and manipulation.

    3. Leverage 3D printing for rapid prototyping and manufacturing, focusing on creating lightweight, modular, and durable components.

Model of the Arm

The robotic arm model used in this project was based on the **DIY Robotics Educative 6-Axis Robot Arm**, which is an educational platform designed to introduce industrial robotics. This model was selected for its versatility and educational value, making it ideal for a project focused on learning robot control and kinematics. 

The robot's mechanical design, including the six degrees of freedom (DOF), is ideal for studying motion planning and robotic kinematics. The arm is actuated using servo motors, and its design allows for easy assembly using 3D-printed components and commonly available hardware.

The complete model, including 3D files for the robot parts and assembly instructions, was sourced from the DIY Robotics community platform, which provides a step-by-step guide to constructing the arm. 

For more information on the original model and instructions, you can visit the [DIY Robotics Educative 6-Axis Robot Arm page]

 

 

Electronics and Control System of the Robot Manipulator

To achieve precise and reliable motion control for the robot manipulator, the electronics design incorporated robust components tailored for the unique requirements of each joint. Here’s an overview of the setup:

Servo Motors

  • Base and Arm Joints (4 DOF) 

    The first four joints, including the base and arm segments, are driven by MG995 servo motors, chosen for their high torque output and stability. These servos are well-suited to handle the load and mechanical stress associated with lifting and positioning the manipulator's arm. 

  • Wrist Joints (2 DOF) 

    The wrist joints, which require precise but less demanding torque, are driven by SG90 micro servos. Their lightweight and compact design make them ideal for these smaller joints. 

Motor Driver and Control

To handle the control of multiple servos simultaneously, a PCA9685 servo driver was integrated into the circuit.

This 16-channel PWM controller allowed precise positioning of all six servos with minimal load on the microcontroller. The key features of the PCA9685 include: 

Microcontroller 

An ESP32 microcontroller serves as the brain of the system.

Its powerful dual-core processor and integrated Wi-Fi capabilities make it an excellent choice for this project

 

 

ROS 2 and MoveIt 2 for the Robotic Arm

To control the robotic arm, we utilize the Robotics Operating System 2nd Version (ROS 2), an open-source framework that supports robot development. Widely used in domains such as autonomous navigation, mapping, and robotic manipulation, ROS 2 facilitates efficient task planning and execution.

For the robotic arm, the MoveIt 2 library serves as the central tool for control and simulation. MoveIt 2 enables seamless integration of inverse kinematics (IK), forward kinematics (FK), motion planning, and path planning, allowing precise manipulation of the arm in three-dimensional environments.

Key Components in ROS 2 Architecture

  1.  
    1.  Robot Description Package:

      This package provides a comprehensive digital representation of the robotic arm, including:

      1. Component Description: Specifications of joints, materials, and physical connections.

      2. 3D Spatial Mapping: A coordinate system for realistic simulations in environments like Gazebo and visualization tools like Rviz.

      3. Coordinate Transformation: Ensures the alignment of digital and physical models.

      4. Command-line Control: Enables efficient joint control through scripting or terminal commands.

    2. MoveIt 2 Integration:

MoveIt 2 orchestrates the robotic arm's movements and ensures task accuracy, encompassing:

  1.  
    1.  
      1. Robot Description File Integration: Imports precise data on the robot's structure.

      2. Motion and Path Planning: Generates optimal trajectories while considering joint constraints and collision avoidance.

      3. Kinematics Solver: Executes FK and IK for precise joint positioning.

      4. Real-world Execution: Translates simulated commands into real-world instructions, ensuring accurate physical operations.

This setup provides a robust framework for developing and testing the robotic arm's capabilities, making it suitable for both simulation and real-world applications.

 

Programming the Robot with MoveIt C++ Interface:

In this section, we will delve into the C++ code snippet provided, explaining the key components and functionalities. The code is responsible for controlling the robotic arm using the Move-It C++ interface, executing a predefined sequence of movements.

#include <rclcpp/rclcpp.hpp>

#include <moveit/move_group_interface/move_group_interface.h>

#include <memory>
 

The code begins by including the necessary libraries, enabling communication with ROS2 and MoveIt.

 void move_to_position(const std::shared_ptr<rclcpp::Node> &node, moveit::planning_interface::MoveGroupInterface &arm_move_group, const std::vector<double> &position)

 

This function, 'move_to_position', is defined to move the robotic arm to a specified joint position. It takes the ROS2 node, the MoveIt 'MoveGroupInterface' for the arm, and the target joint position as parameters.

     bool arm_within_bounds = arm_move_group.setJointValueTarget(position);
 

The function begins by setting the joint values of the robotic arm to the target position. The variable ‘arm_within_bounds’ is a boolean indicating whether the specified joint positions are within the robot's joint limits.

     moveit::planning_interface::MoveGroupInterface::Plan arm_plan;

    bool arm_plan_success = arm_move_group.plan(arm_plan) == moveit::core::MoveItErrorCode::SUCCESS;

A motion planning plan is created, and the `plan()` function is called to compute the trajectory. The variable ‘arm_plan_success’ checks if the planning was successful based on the return value of the planning operation.

     if (arm_plan_success)

    {

        RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Planner Succeed, moving arm and gripper!");

        arm_move_group.move();

        rclcpp::sleep_for(std::chrono::seconds(1)); // Sleep for 1 second

    }

    else

    {

        RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Planner Failed!");

    }

If the planning is successful, it logs a success message, moves the arm using ‘arm_move_group.move()’, and includes a sleep period to ensure stable execution. If planning fails, an error message is logged. 

 void move_robot(const std::shared_ptr<rclcpp::Node> &node)

 

This function, ‘move_robot’, is defined to execute a predefined sequence of movements. It initializes the ‘MoveGroupInterface’ for the robotic arm and specifies several joint positions.

 // Move to pos1

move_to_position(node, arm_move_group, pos1);



// Move to pos2

move_to_position(node, arm_move_group, pos2);



// Move to pos3

move_to_position(node, arm_move_group, pos3);



// Move to pos4

move_to_position(node, arm_move_group, pos4);



// Move to pos5

move_to_position(node, arm_move_group, pos5);



// Move back to home

move_to_position(node, arm_move_group, home);

 

 

The ‘move_robot’ function then calls the ‘move_to_position’ function for each specified joint position, creating a sequence of movements.

 int main(int argc, char **argv)

{

    rclcpp::init(argc, argv);

    std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("simple_moveit_interface");



    move_robot(node);



    rclcpp::spin(node);

    rclcpp::shutdown();

    return 0;

}

 

The “main” function initializes the ROS2 node, calls “move_robot” to execute the predefined movements, enters the ROS2 spin loop, and finally shuts down the node when the program completes.

 

Project Gallery

 

Project information

Flag Counter